(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Building a Map in TurtleBot Simulator

Description: A quick tutorial for how to get SLAM up and running on the TurtleBot in gazebo

Tutorial Level: BEGINNER

Create a Package

Before doing this tutorial you need to install the turtlebot-navigation package, you can do this by entering the following command:

sudo apt-get install ros-<distro>-turtlebot-apps

Replace <distro> with your corresponding ros distribution.

Create a new package and cd into it:

cd ~
mkdir sim_workspace
rosws init ~/sim_workspace /opt/ros/electric
cd ~/sim_workspace
mkdir unversioned
rosws set unversioned --detached
. ~/sim_workspace/setup.bash
cd unversioned
roscreate-pkg turtlebot_gazebo_tutorial turtlebot_gazebo
cd turtlebot_gazebo_tutorial

Next, create a slightly more interesting world file boxes.world with box objects (note that you can lower <updateRate>30</updateRate> to throttle simulation speed to reduce CPU load):

   1 <?xml version="1.0"?>
   2 
   3 <gazebo:world 
   4   xmlns:xi="http://www.w3.org/2001/XInclude"
   5   xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz" 
   6   xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model" 
   7   xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" 
   8   xmlns:window="http://playerstage.sourceforge.net/gazebo/xmlschema/#window" 
   9   xmlns:param="http://playerstage.sourceforge.net/gazebo/xmlschema/#param" 
  10   xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body" 
  11   xmlns:geo="http://willowgarage.com/xmlschema/#geo" 
  12   xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom" 
  13   xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint" 
  14   xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" 
  15   xmlns:ui="http://playerstage.sourceforge.net/gazebo/xmlschema/#ui"
  16   xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering" 
  17   xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable" 
  18   xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
  19   xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics" >
  20 
  21   <thread>4</thread>
  22   <verbosity>5</verbosity>
  23 
  24   <!-- cfm is 1e-5 for single precision -->
  25   <!-- erp is typically .1-.8 -->
  26   <!-- here's the global contact cfm/erp -->
  27   <physics:ode>
  28     <stepTime>0.001</stepTime>
  29     <gravity>0 0 -9.8</gravity>
  30     <cfm>0.0000000001</cfm>
  31     <erp>0.2</erp>
  32     <quickStep>true</quickStep>
  33     <quickStepIters>200</quickStepIters>
  34     <quickStepW>1.0</quickStepW>
  35     <contactMaxCorrectingVel>100.0</contactMaxCorrectingVel>
  36     <contactSurfaceLayer>0.001</contactSurfaceLayer>
  37     <updateRate>300</updateRate> <!-- throttle sim update to 30% real-time -->
  38   </physics:ode>
  39 
  40   <geo:origin>
  41     <lat>37.4270909558</lat><lon>-122.077919338</lon>
  42   </geo:origin>
  43 
  44   <rendering:gui>
  45     <type>fltk</type>
  46     <size>480 320</size>
  47     <pos>0 0</pos>
  48     <frames>
  49       <row height="100%">
  50         <camera width="100%">
  51           <xyz>0.3 0 3</xyz>
  52           <rpy>0 90 90</rpy>
  53         </camera>
  54       </row>
  55     </frames>
  56   </rendering:gui>
  57 
  58 
  59   <rendering:ogre>
  60     <ambient>0.5 0.5 0.5 0.5</ambient>
  61     <sky>
  62       <material>Gazebo/CloudySky</material>
  63     </sky>
  64     <grid>false</grid>
  65     <maxUpdateRate>10.</maxUpdateRate>
  66     <shadowTechnique>none</shadowTechnique>
  67     <shadows>false</shadows>
  68   </rendering:ogre>
  69 
  70   <!-- ground plane -->
  71   <model:physical name="gplane">
  72     <xyz>0 0 0</xyz>    
  73     <rpy>0 0 0</rpy>
  74     <static>true</static>
  75 
  76     <body:plane name="plane">
  77       <geom:plane name="plane">
  78         <laserRetro>2000.0</laserRetro>
  79         <mu1>50.0</mu1>
  80         <mu2>50.0</mu2>
  81         <kp>1000000000.0</kp>
  82         <kd>1.0</kd>
  83         <normal>0 0 1</normal>
  84         <size>51.3 51.3</size>
  85         <segments>10 10</segments>
  86         <uvTile>100 100</uvTile>
  87         <material>Gazebo/GrayGrid</material>
  88       </geom:plane>
  89     </body:plane>
  90   </model:physical>
  91 
  92   <model:physical name="cylinder_1_model">
  93     <xyz>   1.0    0.0    0.0 </xyz>
  94     <rpy>   0.0    0.0   45.0 </rpy>
  95     <body:cylinder name="cylinder_1_body">
  96       <xyz>0 0 0.1</xyz>
  97       <rpy>0 0 0.0</rpy>
  98       <massMatrix>true</massMatrix>
  99       <mass>1.0</mass>
 100       <ixx>0.01</ixx>
 101       <ixy>0.0</ixy>
 102       <ixz>0.0</ixz>
 103       <iyy>0.01</iyy>
 104       <iyz>0.0</iyz>
 105       <izz>0.01</izz>
 106       <cx>0.0</cx>
 107       <cy>0.0</cy>
 108       <cz>0.0</cz>
 109       <geom:cylinder name="cylinder_1_geom">
 110         <xyz>0.0 0.0 0.0</xyz>
 111         <rpy>0.0 0.0 0.0</rpy>
 112         <kp>100000000.0</kp>
 113         <kd>1.0</kd>
 114         <mu1>500.0</mu1>
 115         <mesh>default</mesh>
 116         <size>0.1 0.2</size>
 117         <visual>
 118           <size>0.2 0.2 0.2</size>
 119           <material>Gazebo/LightWood</material>
 120           <mesh>unit_cylinder</mesh>
 121         </visual>
 122       </geom:cylinder>
 123     </body:cylinder>
 124     <static>true</static>
 125   </model:physical>
 126 
 127   <model:physical name="cylinder_2_model">
 128     <xyz>  -0.1   -0.7    0.0 </xyz>
 129     <rpy>   0.0    0.0   45.0 </rpy>
 130     <body:cylinder name="cylinder_2_body">
 131       <xyz>0 0 0.1</xyz>
 132       <rpy>0 0 0.0</rpy>
 133       <massMatrix>true</massMatrix>
 134       <mass>1.0</mass>
 135       <ixx>0.01</ixx>
 136       <ixy>0.0</ixy>
 137       <ixz>0.0</ixz>
 138       <iyy>0.01</iyy>
 139       <iyz>0.0</iyz>
 140       <izz>0.01</izz>
 141       <cx>0.0</cx>
 142       <cy>0.0</cy>
 143       <cz>0.0</cz>
 144       <geom:cylinder name="cylinder_2_geom">
 145         <xyz>0.0 0.0 0.0</xyz>
 146         <rpy>0.0 0.0 0.0</rpy>
 147         <kp>100000000.0</kp>
 148         <kd>1.0</kd>
 149         <mu1>500.0</mu1>
 150         <mesh>default</mesh>
 151         <size>0.1 0.2</size>
 152         <visual>
 153           <size>0.2 0.2 0.2</size>
 154           <material>Gazebo/LightWood</material>
 155           <mesh>unit_cylinder</mesh>
 156         </visual>
 157       </geom:cylinder>
 158     </body:cylinder>
 159     <static>true</static>
 160   </model:physical>
 161 
 162   <model:physical name="box_2_model">
 163     <xyz>  -1.0    0.2    0.0 </xyz>
 164     <rpy>   0.0    0.0    0.0 </rpy>
 165     <body:box name="box_2_body">
 166       <xyz>0 0 0.1</xyz>
 167       <rpy>0 0 0.0</rpy>
 168       <massMatrix>true</massMatrix>
 169       <mass>1.0</mass>
 170       <ixx>0.01</ixx>
 171       <ixy>0.0</ixy>
 172       <ixz>0.0</ixz>
 173       <iyy>0.01</iyy>
 174       <iyz>0.0</iyz>
 175       <izz>0.01</izz>
 176       <cx>0.0</cx>
 177       <cy>0.0</cy>
 178       <cz>0.0</cz>
 179       <geom:box name="box_2_geom">
 180         <xyz>0.0 0.0 0.0</xyz>
 181         <rpy>0.0 0.0 0.0</rpy>
 182         <kp>100000000.0</kp>
 183         <kd>1.0</kd>
 184         <mu1>500.0</mu1>
 185         <mesh>default</mesh>
 186         <size>0.8 0.2 0.2</size>
 187         <visual>
 188           <size>0.8 0.2 0.2</size>
 189           <material>Gazebo/LightWood</material>
 190           <mesh>unit_box</mesh>
 191         </visual>
 192       </geom:box>
 193     </body:box>
 194   </model:physical>
 195 
 196   <model:physical name="box_3_model">
 197     <xyz>   0.2    0.5    0.0 </xyz>
 198     <rpy>   0.0    0.0    0.0 </rpy>
 199     <body:box name="box_3_body">
 200       <xyz>0 0 0.1</xyz>
 201       <rpy>0 0 0.0</rpy>
 202       <massMatrix>true</massMatrix>
 203       <mass>1.0</mass>
 204       <ixx>0.01</ixx>
 205       <ixy>0.0</ixy>
 206       <ixz>0.0</ixz>
 207       <iyy>0.01</iyy>
 208       <iyz>0.0</iyz>
 209       <izz>0.01</izz>
 210       <cx>0.0</cx>
 211       <cy>0.0</cy>
 212       <cz>0.0</cz>
 213       <geom:box name="box_3_geom">
 214         <xyz>0.0 0.0 0.0</xyz>
 215         <rpy>0.0 0.0 0.0</rpy>
 216         <kp>100000000.0</kp>
 217         <kd>1.0</kd>
 218         <mu1>500.0</mu1>
 219         <mesh>default</mesh>
 220         <size>0.9 0.3 0.2</size>
 221         <visual>
 222           <size>0.9 0.3 0.2</size>
 223           <material>Gazebo/LightWood</material>
 224           <mesh>unit_box</mesh>
 225         </visual>
 226       </geom:box>
 227     </body:box>
 228   </model:physical>
 229 
 230   <model:physical name="box_4_model">
 231     <xyz>  -0.8   -0.8    0.0 </xyz>
 232     <rpy>   0.0    0.0  -45.0 </rpy>
 233     <body:box name="box_4_body">
 234       <xyz>0 0 0.1</xyz>
 235       <rpy>0 0 0.0</rpy>
 236       <massMatrix>true</massMatrix>
 237       <mass>1.0</mass>
 238       <ixx>0.01</ixx>
 239       <ixy>0.0</ixy>
 240       <ixz>0.0</ixz>
 241       <iyy>0.01</iyy>
 242       <iyz>0.0</iyz>
 243       <izz>0.01</izz>
 244       <cx>0.0</cx>
 245       <cy>0.0</cy>
 246       <cz>0.0</cz>
 247       <geom:box name="box_4_geom">
 248         <xyz>0.0 0.0 0.0</xyz>
 249         <rpy>0.0 0.0 0.0</rpy>
 250         <kp>100000000.0</kp>
 251         <kd>1.0</kd>
 252         <mu1>500.0</mu1>
 253         <mesh>default</mesh>
 254         <size>0.9 0.3 0.2</size>
 255         <visual>
 256           <size>0.9 0.3 0.2</size>
 257           <material>Gazebo/LightWood</material>
 258           <mesh>unit_box</mesh>
 259         </visual>
 260       </geom:box>
 261     </body:box>
 262   </model:physical>
 263 
 264   <model:physical name="box_5_model">
 265     <xyz>   0.3   -0.8    0.0 </xyz>
 266     <rpy>   0.0    0.0  -20.0 </rpy>
 267     <body:box name="box_5_body">
 268       <xyz>0 0 0.1</xyz>
 269       <rpy>0 0 0.0</rpy>
 270       <massMatrix>true</massMatrix>
 271       <mass>1.0</mass>
 272       <ixx>0.01</ixx>
 273       <ixy>0.0</ixy>
 274       <ixz>0.0</ixz>
 275       <iyy>0.01</iyy>
 276       <iyz>0.0</iyz>
 277       <izz>0.01</izz>
 278       <cx>0.0</cx>
 279       <cy>0.0</cy>
 280       <cz>0.0</cz>
 281       <geom:box name="box_5_geom">
 282         <xyz>0.0 0.0 0.0</xyz>
 283         <rpy>0.0 0.0 0.0</rpy>
 284         <kp>100000000.0</kp>
 285         <kd>1.0</kd>
 286         <mu1>500.0</mu1>
 287         <mesh>default</mesh>
 288         <size>0.1 0.2 0.2</size>
 289         <visual>
 290           <size>0.1 0.2 0.2</size>
 291           <material>Gazebo/LightWood</material>
 292           <mesh>unit_box</mesh>
 293         </visual>
 294       </geom:box>
 295     </body:box>
 296   </model:physical>
 297 
 298 
 299   <!-- White Point light -->
 300   <model:renderable name="point_white">
 301     <xyz>0.0 0.0 8</xyz>
 302     <enableGravity>false</enableGravity>
 303     <light>
 304       <type>point</type>
 305       <diffuseColor>0.5 0.5 0.5</diffuseColor>
 306       <specularColor>.1 .1 .1</specularColor>
 307       <attenuation>0.2 0.1 0</attenuation>
 308       <range>10</range>
 309     </light>
 310   </model:renderable>
 311 
 312 </gazebo:world>

Create robot.launch to bring up default ros nodes for the turtlebot:

   1 <launch>
   2   <param name="robot_description" command="$(find xacro)/xacro.py '$(find turtlebot_description)/urdf/turtlebot.urdf.xacro'" />
   3 
   4   <node name="spawn_turtlebot_model" pkg="gazebo" type="spawn_model" args="$(optenv ROBOT_INITIAL_POSE) -unpause -urdf -param robot_description -model turtlebot" respawn="false" output="screen"/>
   5 
   6   <node pkg="diagnostic_aggregator" type="aggregator_node" name="diagnostic_aggregator" >
   7     <rosparam command="load" file="$(find turtlebot_bringup)/config/diagnostics.yaml" />
   8   </node>
   9   
  10   <node pkg="robot_state_publisher" type="state_publisher" name="robot_state_publisher" output="screen">
  11     <param name="publish_frequency" type="double" value="30.0" />
  12   </node>
  13 
  14 
  15   <!-- The odometry estimator -->
  16 
  17   <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf">
  18     <param name="freq" value="30.0"/>
  19     <param name="sensor_timeout" value="1.0"/>
  20     <param name="publish_tf" value="true"/>
  21     <param name="odom_used" value="true"/>
  22     <param name="imu_used" value="false"/>
  23     <param name="vo_used" value="false"/>
  24     <param name="output_frame" value="odom"/>
  25   </node>
  26 
  27 
  28   <!-- throttling -->
  29   <node pkg="nodelet" type="nodelet" name="pointcloud_throttle" args="load pointcloud_to_laserscan/CloudThrottle openni_manager" respawn="true">
  30     <param name="max_rate" value="20.0"/>
  31     <remap from="cloud_in" to="/camera/depth/points"/>
  32     <remap from="cloud_out" to="cloud_throttled"/>
  33   </node>
  34 
  35   <!-- Fake Laser -->
  36   <node pkg="nodelet" type="nodelet" name="kinect_laser" args="load pointcloud_to_laserscan/CloudToScan openni_manager" respawn="true">
  37     <param name="output_frame_id" value="/camera_depth_frame"/>
  38     <!-- heights are in the (optical?) frame of the kinect -->
  39     <param name="min_height" value="-0.15"/>
  40     <param name="max_height" value="0.15"/>
  41     <remap from="cloud" to="/cloud_throttled"/>
  42   </node>
  43 
  44   <!-- Fake Laser (narrow one, for localization -->
  45   <node pkg="nodelet" type="nodelet" name="kinect_laser_narrow" args="load pointcloud_to_laserscan/CloudToScan openni_manager" respawn="true">
  46     <param name="output_frame_id" value="/camera_depth_frame"/>
  47     <!-- heights are in the (optical?) frame of the kinect -->
  48     <param name="min_height" value="-0.025"/>
  49     <param name="max_height" value="0.025"/>
  50     <remap from="cloud" to="/cloud_throttled"/>
  51     <remap from="scan" to="/narrow_scan"/>
  52   </node>
  53 
  54 
  55 </launch>

Finally, create build_map.launch to start everything needed to build map in simulation:

   1 <launch>
   2   <!-- start gazebo with boxes -->
   3   <param name="/use_sim_time" value="true" />
   4   <node name="gazebo" pkg="gazebo" type="gazebo" args="-u $(find turtlebot_gazebo_tutorial)/boxes.world" respawn="false" output="screen"/>
   5   <include file="$(find turtlebot_gazebo_tutorial)/robot.launch"/>
   6 
   7   <!--- Run gmapping -->
   8   <include file="$(find turtlebot_navigation)/config/gmapping_turtlebot.launch" />
   9 
  10   <!--- Run Move Base  -->
  11   <include file="$(find turtlebot_navigation)/config/move_base_turtlebot.launch" />
  12 
  13 </launch>

Start building a map

To start map building,

roslaunch turtlebot_gazebo_tutorial build_map.launch

You should see turtlebot_boxes.png

See the output

Open a second terminal, setup ROS environment and start rviz with preset mapping views:

. ~/sim_workspace/setup.bash
rosrun rviz rviz -d `rospack find turtlebot_navigation`/nav_rviz.vcg

If you cannot run rviz there are alternative ways to view

Move the robot

In yet another terminal, start the keyboard teleop:

. ~/sim_workspace/setup.bash
roslaunch turtlebot_teleop keyboard_teleop.launch 

After teleoping the turtlebot around a bit, the map should update: turtlebot_map.png

Extensions

Move the TurtleBot using MoveBase

Wiki: turtlebot_simulator/Tutorials/fuerte/Building a Map in TurtleBot Simulator (last edited 2013-08-14 00:11:11 by MarcusLiebhardt)